Skip to content


ai  101  pytorch  classification  nvidia  cuda  install  tensorrt  yolo  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  cmake  gtest  ctest  cpp  c++  format  fmt  multithreading  spdlog  camera  coordinate system  orb  matching  opencv  build  transformation  computer vision  homography  optical flow  of  trackers  cv  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  tips  ign-transport  sensors  lidar  aptly  apt  encryption  pgp  docker  git  bundle  github  hooks  pre-commit  lxd  container  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  snippets  cheat Sheet  python  asyncio  future  click  cli  numpy  project  template  black  isort  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  mock  iterator  generator  logging  tuple  namedtuple  typing  annotation  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  gdb  qos  tag  plugins  msg  node  zero-copy  shm  tutorial  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  rpi  arm  qemu  settings  behavior  plot  visualization  debugging  diagnostic  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  effort  odom  ign  gz  xacro  ros_ign  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  deb  package  setup  local_setup  rosdep  package manager  project settings  vcstool  cross-compiler  nano  texture  tmuxp  rootfs  embedded  zah  linux  rm  ubuntu  ip  ss  network  netstat  snap  deploy  ssh  systemd  mkdocs  extensions  socat  networking  serial  udp  tc  mtu  select  px4  robotics  kalman_filter  kalman  filter  control  todo  vscode-ext  json  yaml  schema  yocto  poky  world  gazebo_ros2_control  position_controller  effort_controller  velocity_controller  urdf  gazebo_ros_force  gazebo_ros_joint_state_publisher  robot_state_publisher  joint_state_publisher  projects  vrx  buoyancy 

ROS2 FastDDS discovery with xml profile


Objective#

  • Show ROS node normal discovery behavior
  • Unicast discovery: Set Node discovery protocol to unicast

For each ROS 2 process running on a computer, one DDS “participant” is created Each DDS participant takes up two unicast ports on the computer.

  • Discovery Unicast port: for discovery / meta-traffic
  • User Unicast port: for user traffic port

ROS2 Node demo#

  • Run Pub/Sub nodes
  • Check open ports
  • Analyze discovery data with wireshark

Domain_ID

Nodes run on domain 0

usage
ros2 run demo_nodes_cpp talker
sudo lsof -i -P -n | grep UDP | grep talker
#
talker    877967            user    9u  IPv4 72699380      0t0  UDP *:7400 
talker    877967            user   10u  IPv4 72699382      0t0  UDP *:7412 
talker    877967            user   12u  IPv4 72699383      0t0  UDP *:7413 
talker    877967            user   14u  IPv4 72699385      0t0  UDP *:60083

The Node/Participant publish multicast discovery data each 3 sec, on port 7400

Multiple node#

terminal1
ros2 run demo_nodes_cpp talker
terminal2
ros2 run demo_nodes_cpp listener

multiple node

if we run more the one node, each of them send multicast discovery data on the the domain port 7400

lsof
sudo lsof -i -P -n | grep UDP | grep 'list\|talker' 
talker    883188            user    9u  IPv4 72872989      0t0  UDP *:7400 
talker    883188            user   10u  IPv4 72872991      0t0  UDP *:7412 
talker    883188            user   12u  IPv4 72872992      0t0  UDP *:7413 
talker    883188            user   14u  IPv4 72872994      0t0  UDP *:34513 
talker    883188            user   15u  IPv4 72872995      0t0  UDP 192.168.1.221:35422 
listener  883200            user    9u  IPv4 72864737      0t0  UDP *:7400 
listener  883200            user   10u  IPv4 72864740      0t0  UDP *:7414 
listener  883200            user   12u  IPv4 72864742      0t0  UDP *:7415 
listener  883200            user   14u  IPv4 72864744      0t0  UDP *:37961 
listener  883200            user   15u  IPv4 72864745      0t0  UDP 192.168.1.221:43254 

Disabled multicast discovery#

To disabled multicast discovery data we need to use fastdds custom profile,
We set the profile by FASTRTPS_DEFAULT_PROFILES_FILE environment variable that point to the profile file

  • The profile disabled multicast discovery
  • Set Node sending discovery unicast data to it’s config peers
usage demo
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/STATIC_profile.xml"
ros2 run demo_nodes_cpp talker

demo#

Run Pub/Talker#

To disabled Node/Participant we need to tale the node where to find the other peer

  • Start nodes on domain_id=0
  • Set the Publisher/Talker node participant number to 20
  • Set the Subscriber/Listener peer node participant number to 22

UNICAST_PROFILE_W.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>20</participantID>
            <builtin>
                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7454</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>
terminal1
source /opt/ros/humble/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/UNICAST_PROFILE_W.xml"
ros2 run demo_nodes_cpp talker
sudo lsof -i -P -n | grep UDP | grep 'list\|talker'
talker    881133            user    9u  IPv4 72808683      0t0  UDP *:7450 
talker    881133            user   10u  IPv4 72808684      0t0  UDP *:7451 
talker    881133            user   12u  IPv4 72808686      0t0  UDP *:56018

We can see that no multicast domain is open, and the node open ports 7450, 7451 according to the domain port calculator

terminal2
source /opt/ros/humble/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/UNICAST_PROFILE_R.xml"
ros2 run demo_nodes_cpp listener

The node send its discovery data to other peer declare at the xml profile in 3 sec interval

for know the peer not running and we got icmp port unreachable message

Running both node#

  • Both node send discovery data in 3 sec interval to each other
sudo lsof -i -P -n | grep UDP | grep 'list\|talker'
talker    881133            user    9u  IPv4 72808683      0t0  UDP *:7450 
talker    881133            user   10u  IPv4 72808684      0t0  UDP *:7451 
talker    881133            user   12u  IPv4 72808686      0t0  UDP *:56018 
talker    881133            user   13u  IPv4 72808687      0t0  UDP 192.168.1.221:42527 
listener  881878            user    9u  IPv4 72822584      0t0  UDP *:7454 
listener  881878            user   10u  IPv4 72822585      0t0  UDP *:7455 
listener  881878            user   12u  IPv4 72822587      0t0  UDP *:51421 
listener  881878            user   13u  IPv4 72822588      0t0  UDP 192.168.1.221:52642 

Profiles#

Publisher/Talker#

UNICAST_PROFILE_W.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>20</participantID>
            <builtin>

                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7454</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>

Subscriber/Listener#

UNICAST_PROFILE_R.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>22</participantID>
            <builtin>
                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7450</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>

Reference#